Note: This tutorial show how to write client for GraspHandleAction action. |
Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags. |
How to write a simple client for opendoors action server
Description: This tutorial shows how to write a simple client for the GraspHandleActionKeywords: move_arm, opendoors, opencupboard
Tutorial Level: INTERMEDIATE
Contents
Code
1 import roslib; roslib.load_manifest('opendoors')
2 import rospy
3 import actionlib
4 import opendoors.msg
5 from geometry_msgs.msg import Pose , PoseStamped
6
7 def main():
8 gripper_client = actionlib.SimpleActionClient('grasp_handle_action',opendoors.msg.GraspHandleAction)
9 print "waiting for server"
10 gripper_client.wait_for_server()
11
12 goal_pose = opendoors.msg.GraspHandleGoal()
13
14 pose_stamped = PoseStamped()
15 pose_stamped.header.frame_id = "torso_lift_link"
16 pose_stamped.header.stamp = rospy.Time.now()
17 pose_stamped.pose.position.x = 0
18 pose_stamped.pose.position.y = 0.7
19 pose_stamped.pose.position.z = 0
20 pose_stamped.pose.orientation.x = 0
21 pose_stamped.pose.orientation.y = 0
22 pose_stamped.pose.orientation.z = 0
23 pose_stamped.pose.orientation.w = 1
24 goal_pose.pose_stamped = pose_stamped
25 goal_pose.arm = "right arm"
26 print "waiting for result"
27 gripper_client.send_goal_and_wait(goal_pose)
28
29 if __name__ == '__main__':
30 rospy.init_node('test_handle_grasp_node')
31 main()
- Now let's break down the code.
These lines are importing things that are necessary for this client.
Here we are creating a node that serves a simple action client for GraspHandleAction and waiting for it to complete initialization.
1 goal_pose = opendoors.msg.GraspHandleGoal()
This is where we create goal which we will subscribe to the action server client we just created. The goal is an GraspHandleGoal and see the specifics at opendoors/GraspHandleGoal.
1 pose_stamped = PoseStamped()
2 pose_stamped.header.frame_id = "torso_lift_link"
3 pose_stamped.header.stamp = rospy.Time.now()
4 pose_stamped.pose.position.x = 0
5 pose_stamped.pose.position.y = 0.7
6 pose_stamped.pose.position.z = 0
7 pose_stamped.pose.orientation.x = 0
8 pose_stamped.pose.orientation.y = 0
9 pose_stamped.pose.orientation.z = 0
10 pose_stamped.pose.orientation.w = 1
11 goal_pose.pose_stamped = pose_stamped
Here we are initializing a PoseStamped for the goal. The position and orientation of the pose was arbitrary but it should be reachable within the frame of reference which was set to "torso_lift_link" in this case. Then we assigns the pose to be a field of the goal we are creating.
1 goal_pose.arm = "right arm"
Here we are setting the goal to take right arm as a field.
1 gripper_client.send_goal_and_wait(goal_pose)
Finally, we are sending the node to the action server client and wait for it for execute the action.